Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Scripting: added VTOL-expo.lua for estimating MOT_THST_EXPO #23701

Open
wants to merge 11 commits into
base: master
Choose a base branch
from

Conversation

tridge
Copy link
Contributor

@tridge tridge commented May 6, 2023

This allows for automatic estimation of MOT_THST_EXPO
Only tested in SITL so far. Expo estimation works well for Callisto model
update: now supports quadplanes as well

libraries/AP_Scripting/applets/VTOL-expo.lua Outdated Show resolved Hide resolved
}

Quaternion q {};
mode_guided.set_angle(q, Vector3f{}, thrust, true);
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I would prefer to add a binding for this full method so it can be used for other things as well.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

the climb_rate_cms_or_thrust is pretty horrible - might be worth trying to come up with a better API

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We can pass const argument in bindings, so we could bind with the true hardcoded and rename to something more useful without having to change copter.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

we could, but I also want bindings that make sense for quadplane. I think we need to think about what guided bindings we want and design a set that are really usable, not just match the current C++ ones for copter, as they are just so weird

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

related to this is the GUID_TIMEOUT hackery, we need a way to set the timeout from scripts properly

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

In general a set_target_attitude_and_thrust() would be more generally useful.

libraries/AP_Scripting/applets/VTOL-expo.lua Outdated Show resolved Hide resolved
@tridge tridge force-pushed the pr-expo-estimator branch 5 times, most recently from bfcd08b to 9b8ec3d Compare May 10, 2023 02:51
@rmackay9
Copy link
Contributor

I've tested this and it's got a small issue with yaw control. The vehicle attempts to face North as it returns to the target location.

@tridge tridge force-pushed the pr-expo-estimator branch 2 times, most recently from 02bbc94 to fa54ba6 Compare May 11, 2023 01:29
if (sitl && is_positive(sitl->vtol_motor_tc.get())) {
const float alpha = calc_lowpass_alpha_dt(1.0 / sitl->loop_rate_hz, 1.0 / sitl->vtol_motor_tc.get());
filtered_command += (command - filtered_command) * alpha;
command = filtered_command;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

We do already slew limit the command up on line 50. Maybe that could be setup to have the desired effect? In any case I think this filtering should be done in the same place as that.

Also we do have the motor test example which allows "virtual" thrust testing, I was planning on using that to match up to real thrust data eventually.

@tridge
Copy link
Contributor Author

tridge commented May 11, 2023

tested on 56kg hybrid hexa from Foxtech:
https://www.youtube.com/watch?v=EHpUuHWWxSU
worked nicely:

2023-05-11 18:27:10.081 Expo: starting tune with expo=0.75
2023-05-11 18:27:17.918 Expo: 0.72 accel=(-2.16,2.47) err=-0.133
2023-05-11 18:27:27.570 Expo: 0.69 accel=(-2.26,2.46) err=-0.095
2023-05-11 18:27:37.850 Expo: 0.67 accel=(-2.13,2.51) err=-0.128
2023-05-11 18:27:47.865 Expo: 0.68 accel=(-2.35,2.64) err=0.040
2023-05-11 18:27:57.716 Expo: 0.68 accel=(-2.25,2.64) err=-0.003
2023-05-11 18:27:57.716 Expo: finished tune 0.68
2023-05-11 18:28:11.882 Expo: saved at 0.68

@tridge tridge force-pushed the pr-expo-estimator branch 2 times, most recently from 3208697 to 2dd56cf Compare May 12, 2023 04:55
this allows simulation of the response time of the VTOL motors to
commands. It appears that real vehicles have response times of the
order of 0.4s
this estimates MOT_THST_EXPO automatically in copter GUIDED mode
when Q_GUIDED_MODE=2 GUIDED mode will start in VTOL if it was in VTOL
when GUIDED is entered. This makes for a much safetr GUIDED mode, so
users don't get fixed wing flight when they don't expect it
get acceleration with no vertical drag
@tridge tridge added DevCallEU and removed WIP labels May 17, 2023
Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

well, I think it's not clear what binding will be best so first one wins.

@tridge tridge removed the DevCallEU label May 17, 2023
@@ -199,8 +199,8 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {

// @Param: GUIDED_MODE
// @DisplayName: Enable VTOL in GUIDED mode
// @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hover at the destination.
// @Values: 0:Disabled,1:Enabled
// @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hhold position while hovering at the destination. If set to 2 then the vehicle will continue hovering if GUIDED mode is entered from a VTOL mode and is hovering. For QRTL and AUTO mode landings it will continue hovering if in the VTOL control part of the landing sequence.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
// @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hhold position while hovering at the destination. If set to 2 then the vehicle will continue hovering if GUIDED mode is entered from a VTOL mode and is hovering. For QRTL and AUTO mode landings it will continue hovering if in the VTOL control part of the landing sequence.
// @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hold position while hovering at the destination. If set to 2 then the vehicle will continue hovering if GUIDED mode is entered from a VTOL mode and is hovering. For QRTL and AUTO mode landings it will continue hovering if in the VTOL control part of the landing sequence.

// @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hover at the destination.
// @Values: 0:Disabled,1:Enabled
// @Description: This enables use of VTOL in guided mode. When enabled the aircraft will switch to VTOL flight when the guided destination is reached and hhold position while hovering at the destination. If set to 2 then the vehicle will continue hovering if GUIDED mode is entered from a VTOL mode and is hovering. For QRTL and AUTO mode landings it will continue hovering if in the VTOL control part of the landing sequence.
// @Values: 0:Disabled,1:Enabled,2:VTOLIfInVTOL
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Maybe "Continue in VTOL"?

@@ -1005,6 +1005,20 @@ void QuadPlane::run_z_controller(void)
last_pidz_init_ms = now;
}
last_pidz_active_ms = now;

#if AP_SCRIPTING_ENABLED
if (thrust_override.start_ms != 0) {
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

If this was above the "last_pidz_active_ms" reset check then you could rely on it to do the reset.

In general I'm not a fan of having this here. The method is called run_z_controller now not only does it not run the Z controller (which we were doing sometimes anyway) it actually runs a different controller. I would prefer to see this in mode_guided.cpp where instead of calling this run_z_controller function it does the throttle override.

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

SITL filter functionality is in the wrong spot (or the existing slew limit is)

I would prefer a new throttle with attitude guided command for more general usefulness.

I would also prefer the new QP functionality to be contained within guided mode.

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

SITL filter functionality is in the wrong spot (or the existing slew limit is)

I would prefer a new throttle with attitude guided command for more general usefulness.

I would also prefer the new QP functionality to be contained within guided mode.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants